Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Contacts - 6D Loop contacts #1309

Open
wants to merge 23 commits into
base: devel
Choose a base branch
from

Conversation

LudovicDeMatteis
Copy link

This PR adds a new type of contact to Crocoddyl.
We defined loop contacts (i.e. between parts of the robot) with 6D constraints (constraint on the contact frames relative position and orientation)

@LudovicDeMatteis LudovicDeMatteis force-pushed the topic/contact-6D-closed-loop branch from cbaace3 to 40327f6 Compare September 24, 2024 15:22
@LudovicDeMatteis LudovicDeMatteis force-pushed the topic/contact-6D-closed-loop branch from 257f608 to 837ac62 Compare October 8, 2024 07:15
@LudovicDeMatteis LudovicDeMatteis force-pushed the topic/contact-6D-closed-loop branch from 837ac62 to edebda5 Compare October 8, 2024 07:16
@@ -399,14 +422,7 @@ void ContactModelMultipleTpl<Scalar>::updateRneaDiff(
assert_pretty(it_m->first == it_d->first,
"it doesn't match the contact name between data and model");
if (m_i->active) {
switch (m_i->contact->get_type()) {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@cmastalli Please have a look here following our discussion

Copy link
Collaborator

@nim65s nim65s left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you provide a test for this, either in C++ or in python ?

@nim65s
Copy link
Collaborator

nim65s commented Oct 8, 2024

An entry in CHANGELOG.md would also be welcome

@LudovicDeMatteis
Copy link
Author

Can you provide a test for this, either in C++ or in python ?

Adding new tests to the factory for these contacts is not direct for me, I will provide a python test for now.

@LudovicDeMatteis
Copy link
Author

I added a Changelog entry, @nim65s let me know if that is enough

Copy link

@Kotochleb Kotochleb left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

calcDiff is still full of memory allocation, being a result of temporary matrices storing the results of multiplications. Those super long operations will have to be split into several smaller ones, but in a somewhat smart way to let compiler properly optimize them. For today, I don't have more time to investigate it and propose some changes, though I will come back to it tomorrow.

For now, it seems ok and seems to be working fine. For the reference, I tested it with Pinocchio v2.7.1.

include/crocoddyl/multibody/contacts/contact-6d-loop.hxx Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/contact-6d-loop.hxx Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/contact-6d-loop.hxx Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/contact-6d-loop.hxx Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/contact-6d-loop.hxx Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/contact-6d-loop.hxx Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/multiple-contacts.hxx Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/multiple-contacts.hxx Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/multiple-contacts.hxx Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/multiple-contacts.hxx Outdated Show resolved Hide resolved
@nim65s
Copy link
Collaborator

nim65s commented Oct 10, 2024

ref. LudovicDeMatteis#2

Copy link

@Kotochleb Kotochleb left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The code looks much better now. The only thing left are dynamic memory allocations

include/crocoddyl/multibody/contacts/contact-6d-loop.hpp Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/contact-6d-loop.hpp Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/contact-6d-loop.hpp Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/contact-6d-loop.hpp Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/contact-6d-loop.hpp Outdated Show resolved Hide resolved
include/crocoddyl/multibody/contacts/contact-6d-loop.hxx Outdated Show resolved Hide resolved
@LudovicDeMatteis
Copy link
Author

@nim65s I added unitests in C++ to the PR. I decided to create a different factory for loop contacts as they are quite different from standard contacts.
I also cherrypicked a commit from Maxime Sabbah's PR to fix an error in updateForce.

@LudovicDeMatteis
Copy link
Author

@Kotochleb most of the code should be fine now, I may have missed or overlook some things though. Let me know if some things should still be changed or if the PR is fine as it is.

@LudovicDeMatteis LudovicDeMatteis force-pushed the topic/contact-6D-closed-loop branch from 4617b2a to 29fbf6e Compare October 11, 2024 22:35
Copy link

@Kotochleb Kotochleb left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Aside from those very minor changes mentioned in this review, everything appears to be all right. I ran unittests for the code compiled in both Release with -O3 and Release with -O3 -march=native -mavx -mfma. Both cases are passing. The same goes for dynamic memory allocation and and matrix resizing checks from Eigen. If the suggestions will be resolved I will approve the PR

Remove bindings for old data and change operation order for dvel_dq
@LudovicDeMatteis
Copy link
Author

Aside from those very minor changes mentioned in this review, everything appears to be all right. I ran unittests for the code compiled in both Release with -O3 and Release with -O3 -march=native -mavx -mfma. Both cases are passing. The same goes for dynamic memory allocation and and matrix resizing checks from Eigen. If the suggestions will be resolved I will approve the PR

I made these changes @Kotochleb. I compiled in Debug just fine

@cmastalli cmastalli assigned cmastalli and unassigned cmastalli Nov 5, 2024
@cmastalli cmastalli self-requested a review November 5, 2024 10:17
Copy link
Member

@cmastalli cmastalli left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

First of all, thanks for pushing this relevant feature, @LudovicDeMatteis!

This PR handles closed-loop kinematics based on an implicit method, which certainly looks like our acceleration-based scleronomic contact constraints. However, there are small, yet important differences, i.e.,

  • "Closed-loop kinematics (or a chord) produces constraint forces in two bodies"

Moreover, in a general connectivity graph, we have a cluster composed of more than one close-loop kinematics (or chords). Each chord can be defined by two bodies that are constrained, with forces that, of course, propagate in each of them.

In short, I propose extending these notions to our "contact abstract class". To simplify the changes, I describe the action task for the simple case of a cluster with a single chord (your work) below. But, perhaps, we should later make it better. Let's discuss this in a meeting.

  1. Rename ContactModelAbstractTpl to KinematicConstraintModelAbstractTpl and ContactDataAbstractTpl to KinematicConstraintDataAbstractTpl. This involves a deprecation procedure for the ContactModelAbstractTpl and ContactDataAbstractTpl.
  2. Rename ContactItemTpl to KinematicConstraintItemTpl. This includes the deprecation of ContactItemTpl.
  3. Rename ContactModelMultipleTpl to KinematicConstraintModelMultipleTpl and ContactDataMultipleTpltoKinematicConstraintDataMultipleTpl. Again, it involves a deprecation procedure for ContactModelMultipleTplandContactDataMultipleTpl`
  4. Update unit test given changes in 1, 2, 3, and 4. This includes renaming files.
  5. Introduce a std::list for the two bodies' frame IDs and placements in https://github.com/loco-3d/crocoddyl/blob/devel/include/crocoddyl/multibody/contact-base.hpp#L174-L175. This involves adapting setter and getter functions. Note that it assumes a single chord per cluster.
  6. Introduce the notion of a list of forces in ForceDataAbstractTpl. This will allow us to store fext for the two bodies. To do this, our KinematicConstraintModelAbstract needs to include the notion of "the number of constrained forces".
  7. Introduce a std::list for a0 and da0_dx for each body in https://github.com/loco-3d/crocoddyl/blob/devel/include/crocoddyl/multibody/contact-base.hpp#L212-L213. Optionally, we could take the opportunity to rename a0 and da0_dx to ac and dac_dx, respectively.
  8. Rename ContactModel6DLoopTpl to KinematicLoopModelTpl. Same for the data structure.
  9. Simplify ContactModel6DLoopTpl and ContactData6DLoopTpl by reusing the objects in the KinematicConstraintModelAbstractTpl, ForceDataAbstractTpl, and KinematicConstraintDataAbstractTpl classes. This requires changes in the Python bindings.

Unfortunately, I am asking for a bunch of painful things to develop. I am sorry about this and am open to discussing possibilities. However, I must say that this type of work should be done together to avoid these types of "extreme" changes.

I thank you for your effort, @LudovicDeMatteis and @nmansard! I am really interested in having such a feature in Crocoddyl, as you guys do. But, I believe we need to do it better.

I'll be in humanoids, perhaps we can also further discussing this topic there

ContactModel6DLoopTpl(boost::shared_ptr<StateMultibody> state,
const int joint1_id, const SE3 &joint1_placement,
const int joint2_id, const SE3 &joint2_placement,
const pinocchio::ReferenceFrame ref,
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

To be consistent with other contacts, let's rename this to type, e.g.,

Suggested change
const pinocchio::ReferenceFrame ref,
const pinocchio::ReferenceFrame type,

Please adapt the documentation, other constructors, and Python bindings appropriately.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Keeping this for the discussion for now

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Following last week discussion, I changed ref to type to remain consistent with other contacts API. If we need some renaming, this should be done in another PR for refactoring

Comment on lines 65 to 76
pinocchio::updateFramePlacements<Scalar>(*state_->get_pinocchio().get(),
*d->pinocchio);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is very inefficient. We should update the frame placements for joints 1 and 2.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I removed this since we actually didn't need frame placements (but only joint placements)

Comment on lines 67 to 78
d->j1Xf1.noalias() = joint1_placement_.toActionMatrix();
d->j2Xf2.noalias() = joint2_placement_.toActionMatrix();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We are not interested in storing these values, but their inverses. Moreover, their inverses are constant and should be computed when creating data. See this example: https://github.com/loco-3d/crocoddyl/blob/devel/include/crocoddyl/multibody/contact-base.hpp#L193

As a final note, we are not using id or fXj from the base class. We should pick the joint 1 to store these values, similar spirit to the development in the paper. This indeed leads to many other comments such as

  • We should use get/set_reference and get/set_id to store joint 1 information.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Indeed, I changed the way values are stored and computed. For the final note, I suggest that we wait for the discussion in case anything changes on that.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Adding a comment for the final note. As discussed, we are using parent joint id and relative placement to identify the contact points here. However, Base::id is a FrameIndex not a jointIndex, so it cannot be used directly. I suggest we wait for a larger refactoring to change this properly.

gains_[1] *
(joint1_placement_.toActionMatrixInverse() * d->v1_partial_dq -
d->f1Mf2.act(d->f2vf2).toActionMatrix() *
(d->f1Jf1 - d->f1Xf2 * d->f2Jf2) -
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is inefficient. We should use Jc.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This comment is on outdated code, it has been changed since

d->f1Xf2 * joint2_placement_.toActionMatrixInverse() *
d->v2_partial_dq);
d->da0_dx.rightCols(nv).noalias() +=
gains_[1] * (d->f1Jf1 - d->f1Xf2 * d->f2Jf2);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same here, let's use Jc.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same here, the code is outdated

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants